Skip to content


tag  jupyter  tips  ai  deep learning  beginner  regression  reinforcement learning  q learning  gym  gymnasium  ardupilot  None  ros2  dds  micro ros  xrce  sitl  plugin  SITL  debug  rangefinder  pymavlink  mavros  gazebo  distance sensor  system_time  timesync  garden  cmake  gtest  ctest  101  cpp  c++  format  fmt  multithreading  spdlog  cyclonedds  eprosima  fastdds  simulation  config  ignition  bridge  sdf  ign-transport  camera  sensors  lidar  aptly  apt  repository  repo  local  mirror  encryption  pgp  docker  container  state  networking  network  nvidia  python  app  devcontainer  gui  tutorial  volume  mount  compose  multi-stage  stage  docker compose  git  bundle  submodules  github  hooks  pre-commit  lxd  lxc  x11  profile  vscode  marpit  presentation  marp  markdown  mermaid  mkdocs  video  ffmpeg  gstreamer  cheat-sheet  sdp  v4l2loopback  gi  kml  geo  gis  spatial  gdal  ogr  raster  vector  snippets  cheat Sheet  asyncio  future  click  cli  cupy  numpy  gpu  dev container  deb  debian  package  setup  stdeb  project  hydra  yaml  configuration  matplotlib  3d  subplot  template  black  isort  templates  cookiecutter  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  from a-z  fixture  scope  logging  pytest.ini  mock  enum  flag  iterator  generator  yml  logging config  tuple  namedtuple  typing  annotation  generic  literal  protocol  self  typed dict  typevar  pyzmq  zmq  msgpack  action  namespace  remap  control2  ros2_control  effort  velocity  gdb  qos  plugins  msg  node  zero-copy  shm  algorithm  calibration  diff  pid  dev  colcon  colcon_cd  settings  behavior  py_trees  bt  behavior_trees  blackboard  plot  visualization  debugging  diagnostic  DiagnosticTask  diagnostics  tutorials  gst  math  apm  rat_runtime_monitor  bag  rosbag  rosbags  tools  ros  web  rosbridge  vue  binding  discovery  gazebo-classic  launch  spawn  model  cook  gps  imu  ray  gazebo_ros_ray_sensor  ultrsonic  range  ultrasonic  gazebo classic  wrench  odom  gz  world  vscode tips  ign  xacro  diff_drive  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  nav  slam  test  rclpy  goal abort  cancel goal  action client  action server  custom messages  executor  MultiThreadedExecutor  SingleThreadedExecutor  param  dynamic-reconfigure  service  client  setup.py  package.xml  parameter  parameters  custom  msgs  executers  pub  sub  rqt  rviz  rviz2  pose  marker  tf2  local_setup  rosdep  package manager  project settings  vcstool  urdf  robot_state_publisher  urdf_to_graphiz  joint  link  zenoh  tags  hands on  webinar  cross-compiler  nano  rpi  texture  joints  tmuxp  loop device  rootfs  embedded  zah  linux  rm  ubuntu  sudo  sudoers  nopasswd  visudo  udev  key  gpg  sign  commands  update-alternative  dpkg  ip  ss  netstat  snap  deploy  ssh  systemd  socat  serial  udp  tc  mtu  select  robotics  path planning  trajectory  speed  kalman_filter  kalman  filter  control  code  extensions  json  schema  yocto  poky  qemu  projects  courses to follow  matrix  graphics  rotation  2d  drone  quad  uav  design  vrx  buoyancy 

Table of Content

ros2_shm_demo/
├── CMakeLists.txt
├── LICENSE
├── msg
│   └── ShmTopic.msg
├── package.xml
└── src
    ├── listener.cpp
    └── talker.cpp

msg#

ShmTopic.msg
# A generic char array allows passing arbitrary data.
#
char[256] data
uint8 size
uint64 counter

uint8 MAX_SIZE=255

src#

talker#

talker.cpp
#include <chrono>
#include <cstring>
#include <memory>
#include <string>
#include <utility>

#include "rclcpp/rclcpp.hpp"

#include "ros2_shm_demo/msg/shm_topic.hpp"

using namespace std::chrono_literals;

class Talker : public rclcpp::Node {
private:
  using Topic = ros2_shm_demo::msg::ShmTopic;

public:
  explicit Talker(const rclcpp::NodeOptions &options)
      : Node("shm_demo_talker", options) {

    auto publishMessage = [this]() -> void {
      auto loanedMsg = m_publisher->borrow_loaned_message();

      populateLoanedMessage(loanedMsg);

      m_publisher->publish(std::move(loanedMsg));
      m_count++;
    };

    rclcpp::QoS qos(rclcpp::KeepLast(10));
    m_publisher = this->create_publisher<Topic>("chatter", qos);
    m_timer = this->create_wall_timer(1s, publishMessage);
  }

private:
  uint64_t m_count = 1;
  rclcpp::Publisher<Topic>::SharedPtr m_publisher;
  rclcpp::TimerBase::SharedPtr m_timer;

  void populateLoanedMessage(rclcpp::LoanedMessage<Topic> &loanedMsg) {
    Topic &msg = loanedMsg.get();

    // Create the data.
    // In general this will not be constant.
    // Ideally we would create it in place but the ROS API does not allow
    // that. Therefore we need to copy it to the loaned message.

    std::string payload{"Hello World"};

    // We can track a quasi dynamic (bounded) size like this to avoid
    // copying more data than needed.
    msg.size = (uint8_t)std::min(payload.size(), (size_t)Topic::MAX_SIZE);
    msg.counter = m_count;

    // Note that msg.data is a std::array generated by the IDL compiler
    std::memcpy(msg.data.data(), payload.data(), msg.size);

    RCLCPP_INFO(this->get_logger(), "Publishing %s %lu", payload.c_str(),
                msg.counter);
  }
};

int main(int argc, char *argv[]) {
  rclcpp::init(argc, argv);
  rclcpp::NodeOptions options;
  rclcpp::spin(std::make_shared<Talker>(options));
  rclcpp::shutdown();

  return 0;
}

listener#

listener.cpp
#include <cstring>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "ros2_shm_demo/msg/shm_topic.hpp"

class Listener : public rclcpp::Node {
private:
  using Topic = ros2_shm_demo::msg::ShmTopic;

public:
  explicit Listener(const rclcpp::NodeOptions &options)
      : Node("shm_demo_listener", options) {

    // subscription callback to process arriving data
    auto callback = [this](const Topic::SharedPtr msg) -> void {
      // Read the message and perform operations accordingly.
      // Here we copy the data and display it.

      std::memcpy(m_lastData, msg->data.data(), msg->size);
      m_lastData[Topic::MAX_SIZE] =
          '\0'; // in case there was no zero termination

      RCLCPP_INFO(this->get_logger(), "Received %s %lu", m_lastData,
                  msg->counter);
    };

    rclcpp::QoS qos(rclcpp::KeepLast(10));
    m_subscription = create_subscription<Topic>("chatter", qos, callback);
  }

private:
  rclcpp::Subscription<Topic>::SharedPtr m_subscription;

  char m_lastData[256];
};

int main(int argc, char *argv[]) {
  rclcpp::init(argc, argv);
  rclcpp::NodeOptions options;
  rclcpp::spin(std::make_shared<Listener>(options));
  rclcpp::shutdown();

  return 0;
}

CMakeLists#

cmake_minimum_required(VERSION 3.8)
project(ros2_shm_demo)
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(rclcpp REQUIRED)

include_directories(include)
#msg
set(msg_files
  "msg/ShmTopic.msg"
)

rosidl_generate_interfaces(${PROJECT_NAME}
  ${msg_files}
)
ament_export_dependencies(rosidl_default_runtime)

# talker
add_executable(talker
   src/talker.cpp
)
ament_target_dependencies(talker
   "rclcpp"
)
rosidl_get_typesupport_target(cpp_typesupport_target "${PROJECT_NAME}" "rosidl_typesupport_cpp")
target_link_libraries(talker
  ${cpp_typesupport_target}
)
install(TARGETS talker DESTINATION lib/${PROJECT_NAME})

# listener
add_executable(listener
  src/listener.cpp
)

ament_target_dependencies(listener
  "rclcpp"
)
rosidl_get_typesupport_target(cpp_typesupport_target "${PROJECT_NAME}" "rosidl_typesupport_cpp")
target_link_libraries(listener
  ${cpp_typesupport_target}
)
install(TARGETS listener DESTINATION lib/${PROJECT_NAME})

endif()

ament_package()